-
Notifications
You must be signed in to change notification settings - Fork 17.9k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
AP_ExternalControl: initial implementation of external control library #24549
Conversation
4d61d20
to
c6a18da
Compare
/* | ||
set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw | ||
velocity is in earth frame, NED, m/s | ||
*/ |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Should also say the frame convention for yaw rate? Even @lthall has realized the mavlink API's are not quite cut and dry. Although I don't recommend reading too much of this thread, this comment is useful.
mavlink/mavlink#2013 (comment)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Yeh, I am going to put a PR in to fix this mistake. Once I saw it I wonder why I missed it the first time.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Nice. Please tag me, so we can follow the same convention here.
libraries/AP_DDS/AP_DDS_Client.cpp
Outdated
Vector3f linear_velocity { | ||
float(rx_velocity_control_topic.twist.linear.y), | ||
float(rx_velocity_control_topic.twist.linear.x), | ||
float(-rx_velocity_control_topic.twist.linear.z) }; | ||
const float yaw_rate = -rx_velocity_control_topic.twist.angular.z; | ||
external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Here are the test results for the frame orientations:
Positive x (correctly went East):
Positive y (correnctly went North):
Negative z (Wrongfully went Up):
Positive Yaw (correctly went CounterClockwise looking from above):
Thus, simply changing the linear z axis should solve it.
Vector3f linear_velocity { | |
float(rx_velocity_control_topic.twist.linear.y), | |
float(rx_velocity_control_topic.twist.linear.x), | |
float(-rx_velocity_control_topic.twist.linear.z) }; | |
const float yaw_rate = -rx_velocity_control_topic.twist.angular.z; | |
external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate); | |
Vector3f linear_velocity { | |
float(rx_velocity_control_topic.twist.linear.y), | |
float(rx_velocity_control_topic.twist.linear.x), | |
float(rx_velocity_control_topic.twist.linear.z) }; | |
const float yaw_rate = -rx_velocity_control_topic.twist.angular.z; | |
external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Also tested to see if the frame orientations were consistent with #23541. Everything except the z linear axis is perfect
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Here are the test results for the frame orientations: Positive x (correctly went East): Positive y (correnctly went North): Negative z (Wrongfully went Up): Positive Yaw (correctly went CounterClockwise looking from above):
Thus, simply changing the linear z axis should solve it.
This negative for Z should go in the copter API. The external AHRS said positive Z is down, and copter implements it differently.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This negative for Z should go in the copter API. The external AHRS said positive Z is down, and copter implements it differently.
Yes, we should definatly be using NED where positive Z is down. It can get a bit mixed up because positive altitude is up and I have not converted the position controller to NED yet but I have done most of the work in the background to make that happen. I intend it to be done by the time we fix the units.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The suggestion from Pedro would solve it for Copter but break other vehicles. I have added a negative in the Copter implementation in this commit, as well as a comment why.
b4251a1
If/When copter transitions to NED for velocity control, the interface in AP_ExternalControl will not change, because it's already NED.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@pedro-fuoco In my testing, I see positive X going west.
c6a18da
to
657d9da
Compare
After taking a deeper review:
|
bc92988
to
8185ba6
Compare
After some discussion with @lthall and Steve (lead of ROS2 navigation framework), and reading REP147, we're put in an interesting position.
Given these conflicts, we decided the following is a best approach for the first PR:
|
} | ||
|
||
|
||
#endif // AP_DDS_ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Missing newline.
7d4f687
to
f5f491b
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Just re-tested everything with the ros2 cli. ENU is being followed perfectly and it is nice to filter the messages by frame_id (in this case, ignoring everything that isn't "map" frame). It will make the body-frame version of this easier to implement.
The command I used to test it was:
ros2 topic pub /ap/cmd_vel geometry_msgs/msg/TwistStamped '{header: {frame_id: "map"}, twist: {linear: {x: 1}}}'
LGTM!
ac46597
to
d5b1ef9
Compare
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com> Co-authored-by: Andrew Tridgell <tridge60@gmail.com>
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com> Co-authored-by: Andrew Tridgell <tridge60@gmail.com>
d5b1ef9
to
38a796d
Compare
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com> Co-authored-by: Andrew Tridgell <tridge60@gmail.com>
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
38a796d
to
b9afe37
Compare
This is a very basic implementation of an external control library, just to unblock @pedro-fuoco
Relates to #23363
Testing Instructions
Run sim_vehicle with --enable-dds --console --map
Set DDS_ENABLED param to 1
Use mavproxy to arm the vehicle, set the mode to guided, and takeoff to ~50m
Run the microROS agent like normal
Verify with ros2 CLI that you see the
ap/cmd_vel
topicPublish commands to
ap/cmd_vel
, or use rqt. Current behavior is thisWe do need to decide if the cmd_vel topic should be in body frame or map frame. According to REP-147, the cmd_vel topic i in body frame. Perhaps we should use the frame ID to either
body
ormap
for these different ones? Or a different topic? We have to decide based on clarity (topics are easier to notice than frame ID's), but additional subscribers impact flash, code size, and RAM/CPU usage. https://ros.org/reps/rep-0147.html#rate-interface